(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Sharing Resources Between Different State Editors

Description: Shows you how to share system resources between different state editors through run_rcommander's robot parameter.

Tutorial Level: INTERMEDIATE

Next Tutorial: Simplifying Integration of ROS Actions with SimpleStateBase

Why share resources between different state editors?

In this mini-tutorial, we will discuss sharing resources between different State editors in RCommander. Frequently in ROS we will need to initialize various network clients to communicate to other parts of our system and it would be more efficient, or even necessary, to share those resources rather than reinitializing them in each state editor. RCommander facilitates this by taking in a generic object instance and will pass it to any state that declares a set_robot method.

Creating a Shared Object

We begin by modifying our standard RCommander initialization file from the previous tutorials (my_rcommander.py):

   1 import roslib; roslib.load_manifest('my_rcommander')
   2 import rcommander.rcommander as rc
   3 import rospy
   4 import tf
   5 
   6 class MyRobotClass:
   7     def __init__(self):
   8         self.some_resource = "hello"
   9 
  10 rospy.init_node('my_rcommander', anonymous=True)
  11 robot = MyRobotClass()
  12 rc.run_rcommander(['default', 'myrobot'], robot)

Here, the change from the basic initialization is the addition of a robot parameter to the run_rcommander method. To use this new resource in our states open my_sleep_tool.py and insert the set_robot method below into MySleepSmachState.

   1 import smach
   2 import rospy
   3 
   4 class MySleepSmachState(smach.State):
   5 
   6     def __init__(self, sleep_time):
   7         smach.State.__init__(self, outcomes=['preempted', 'done'], input_keys=[], output_keys=[])
   8         self.sleep_time = sleep_time
   9 
  10     def execute(self, user data):
  11         #Use our new resource!
  12         print 'Using', self.robot.some_resource, '!'
  13         r = rospy.Rate(30)
  14         start_time = rospy.get_time()
  15         while (rospy.get_time() - start_time) < self.sleep_time:
  16             r.sleep()
  17             if self.preempt_requested():
  18                 self.services_preempt()
  19                 return 'preempted'
  20         return 'done'
  21 
  22     def set_robot(self, robot):
  23         self.robot = robot

In the above, robot is just simply the object that we passed to run_rcommander. You now have the basics of creating new capabilities in RCommander, congratulations! However, if you want to be a TRUE expert, proceed to the next tutorial: Simplifying Integration of ROS Actions with SimpleStateBase.

Wiki: rcommander_core/tutorials/Sharing Resources Between Different States Editors (last edited 2012-04-16 16:49:57 by HaiDNguyen)